Collision Meshes for simulating robots in Gazebo

Adam Conkey
7 min readJan 16, 2021

This is a step-by-step guide for processing mesh files in MeshLab for real-time simulation in Gazebo. You can find all meshes, URDFs, and associated files in my GitHub repo.

The Problem

Most mesh resources you can get your hands on (e.g. generated from CAD models, 3D Warehouse, etc.) look nice, but are problematic for physics simulators. The models often include intricate features and complex geometries that are a nightmare for modeling contact dynamics. Let’s look at the KUKA iiwa robot in Gazebo:

KUKA iiwa in Gazebo using visual meshes as collision meshes (real-time factor is 0.02)

Here I am using the same visual models that you see as the collision models. Take note of the real-time factor highlighted in yellow. The real-time factor tells you how fast the simulation is stepping in time relative to how things would behave in the real world. A value of 1.0 means the simulation is running just like you would experience it in the real world, a value in the range [0.0, 1.0) means it is running slower than real-time, and a value greater than 1.0 means it is in super-realtime. Using the visual meshes as collision models, we are at 0.02. That, is abysmal. We can do better.

Preliminaries

If you want to run this on your own machine, you’ll need to make sure a few things are installed first. If you’re just reading the text and looking at the pretty pictures, feel free to skip ahead to the next section.

I’m going to assume you have some basic familiarity with ROS and building catkin workspaces. I also assume you’re on Ubuntu 18.04 and ROS Melodic. Here are some apt installs:

sudo apt install meshlab ros-melodic-desktop ros-melodic-gazebo11-ros ros-melodic-gazebo11-ros-control

Note that Gazebo11 is important if you want to use the DART physics engine, which I strongly recommend. The contact dynamics for manipulation are much, much better in DART than the ODE default. DART comes included in Gazebo11 now so you don’t have to build from source.

You can then clone the GitHub repo into a catkin workspace (the following assumes it’s called catkin_ws and located in your home directory) and build it:

cd $HOME/catkin_ws/src
git clone https://github.com/adamconkey/blog.git
catkin build
source $HOME/catkin_ws/devel/setup.bash

All of the relevant files are in blog/robots_description.

Making Better Collision Models

We’ll use MeshLab to edit the meshes. There are likely better mesh editing programs, but I’ve come to rely on MeshLab because it’s free, works well on Ubuntu, and performs every operation I’ve ever needed to do. Let’s look first at the base link of the robot:

roscd robots_description/meshes/iiwa/visual
meshlab link_0.stl
Original visual mesh for the base link of the KUKA iiwa robot in MeshLab

If you look at the bottom of the base link, you’ll see the mount points for the robot are raised and the features are relatively detailed:

Bottom view of base link in MeshLab

While it is accurate from a modeling perspective, it is bad for simulation! Let’s look at the contacts rendered in Gazebo.

roslaunch robots_description bad_iiwa.launch
Contacts of base link rendered in Gazebo

Each blue ball is a contact, and the green lines show the force vector active at each contact. The detailed features in the mesh around the mount points are causing an unusual number of contacts being rendered. This is the primary reason why the real-time simulation factor has tanked to a near standstill. This is particularly silly, because it’s a fixed joint between the robot and the world — it’s never going to move from that spot! Let’s fix it.

The first thing we’ll do is take the convex hull of the mesh. This will get rid of all the intricacies of the mesh complicating the contact dynamics. In MeshLab, select Filters > Remeshing, Simplification and Reconstruction > Convex Hull. We get the following:

Convex hull of base link from top view (left) and bottom view (right)

To save the mesh, select File > Export Mesh As… and select the path. In my case this is robots_description/meshes/iiwa/collision/link_0.stl. If we look at the contacts in Gazebo again, we can see things have improved:

Gazebo contacts using convex hull for collision model of base link

Note there are far fewer contacts than before, and the real-time factor has gone up to 0.71. Pretty good! But, we can do even better.

If you look at the bottom panel in MeshLab, it tells you how many faces the mesh has. The convex hull mesh at this point has 716 faces. That’s not unreasonable, and a great improvement over the nearly 10,000 faces it had originally, but for such a simple geometry it’s still excessive. We can reduce the number of faces by selecting Filters > Remeshing, Simplification and Reconstruction > Simplification: Quadratic Edge Collapse Decimation. This will bring up a popup like this:

As a guiding principle, you want to set Target number of faces as low as you can while still maintaining the geometry of the object. I usually find 100 to be a good target to try, though for this link you could likely get away with fewer. Once you set the target number of faces, click Apply and then Close. The mesh with 100 faces looks like this:

Base link mesh with 100 faces

You can see it still retains the basic geometry of the link but now has 100 faces, compared to the nearly 10,000 faces our original visual mesh had. The real question is, did it help our simulation? Well:

Gazebo contacts for base link using simplified collision model

You can see the number of contacts has reduced dramatically, AND, check out that real-time factor. We’re at 1.0! With just a couple mesh manipulations we went from watching paint dry to a real-time simulation.

We only modified the base link mesh so far, but similar issues will arise with the other links as soon as they come in contact with something in the environment. A similar procedure can be used for the remaining links, giving the following results:

Visual and collision meshes for all links
Full collision model in rviz

It’s not as attractive as using the visual meshes, but simulating collision dynamics with this model is far easier, and the end result is a much faster simulation in Gazebo. And they don’t need to be pretty! You will only see the visual models in the visual simulation rendering while the collision models are used for the backend contact modeling.

Extra Tips

Sometimes you can get some weird artifacts when doing face reduction:

Face reduction artifact

If that happens, I’ve found two helpful things. First, you can flip the order of operations and first do a face reduction, then convex hull. You may end up with a mesh that doesn’t fully encapsulate the visual model if your face reduction is aggressive, but you’ll end up with something close. I had to do this flipped procedure for some of the intermediate meshes. Another trick is to do one extra simplification step before face reduction. Select Filters > Remeshing, Simplification and Reconstruction > Simplification: Clustering Decimation. You should see a window like this:

I just took the default options and hit Apply and then Close. This results in a smoother mesh like this:

Mesh after clustering decimation

Now the face reduction procedure can be applied and hopefully the strange artifacts are gone.

There are likely some other helpful operations in MeshLab. If you’re struggling to get a nice collision mesh, it may be worth just trying different operations with their default values and see what the outcome is (that is, after all, how I figured out the procedure I described). One unfortunate thing about MeshLab is there doesn’t seem to be an undo feature! When I make a mistake or don’t like the outcome, I just exit out and start over without saving the mesh.

Final Thoughts

I used both convex hull and face reduction in part to show the impact of each. Convex hull can help the simulation somewhat, as we saw with the base link, but in the end the number of faces will have a great impact. You could skip the convex hull step altogether and end up with some nice collision models, or maybe you just take the convex hull. It all depends on the complexity and quality of your initial model.

The collision models we ended up with are suitable for a robot arm because in many robotics applications it’s desirable to avoid collisions. That means we are unlikely to be performing many dexterous manipulations with the arm itself, and we can get away with a somewhat boxy over-conservative collision model. However, if you are processing collision models for an end-effector like a gripper or multi-fingered hand, you want to ensure your mesh simplification stays true to the original mesh geometry so manipulations behave as you expect. The same is true for processing objects in the environment that you want to manipulate. There is a balance to strike between collision models with really simple contact dynamics for fast simulation, and sufficiently complex models that allow realistic interactions.

--

--

Adam Conkey

PhD student interested in robotics, AI, machine learning, and reinforcement learning. adamconkey.github.io